Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add new joint range limiter for hardware interfaces #5

Open
wants to merge 41 commits into
base: add-simple-joint-limiter
Choose a base branch
from

Conversation

saikishor
Copy link

Add new hardware joint range limiter to integrate in the resource_manager

Copy link

@destogl destogl left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I was going the same way with JointStaturation Limiter when extending for double limits. What I see here that we have very similar calculation in the RangeLimmiter and the JointSaturationLimiters. So here the question. Why not to add additional on_enfoce method to the interface that implements also this kind of limiting and then extend JointSatutrationLimiter (where we reuse most of the calculations).

This way we make sure that when we implement actually another type of limiter, we will make sure that all methods are implemtend too.

@@ -70,55 +69,58 @@ class JointLimiterInterface
// TODO(destogl): get limits from URDF

// Initialize and get joint limits from parameter server
for (size_t i = 0; i < number_of_joints_; ++i)
if (has_parameter_interface())
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why to check this? is it possible that this happens? This is a mandatory paramter, so I would propose to check this differently, i.e., not add big if, but just exit the method with error if this argument is not correct.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we are integrating this inside the ResourceManager/ResourceStorage right now we don't have this, and may be we don't want to log things in realtime, that's one more reason for it to check if this interface is set or not. I think it is important.

node_logging_itf_ = logging_itf;
updated_limits_.writeFromNonRT(joint_limits_);

if ((number_of_joints_ != joint_limits_.size()) && has_logging_interface())
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we should check if logger is provided differently. This is a bit strange way to do that. Maybe to add setter that returns error if value is not correct. Because we are checking function arguments using external method. I don't find this very nicely solved.

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

And also you are doing check after everyting is assigned. Should't we do this at the begin of the method?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I can change it to use it properly. This is a new init method and this will take a vector of LimitsType and you will need to check if this size is good or not w.r.t joint_names size

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's add the JointLimits into the SoftLimits

* \param[in,out] desired_joint_states physical quantity that should be adjusted to obey the
* limits. \returns true if limits are enforced, otherwise false.
*/
JOINT_LIMITS_PUBLIC bool on_enforce(std::vector<double> & /*desired_joint_states*/) override;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

here we shouldn't have the argument name commented out.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK make sense. I will remove it

Copy link

@destogl destogl left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I was going the same way with JointStaturation Limiter when extending for double limits. What I see here that we have very similar calculation in the RangeLimmiter and the JointSaturationLimiters. So here the question. Why not to add additional on_enfoce method to the interface that implements also this kind of limiting and then extend JointSatutrationLimiter (where we reuse most of the calculations).

This way we make sure that when we implement actually another type of limiter, we will make sure that all methods are implemented too.

@saikishor
Copy link
Author

saikishor commented Apr 10, 2024

I was going the same way with JointStaturation Limiter when extending for double limits. What I see here that we have very similar calculation in the RangeLimmiter and the JointSaturationLimiters. So here the question. Why not to add additional on_enfoce method to the interface that implements also this kind of limiting and then extend JointSatutrationLimiter (where we reuse most of the calculations).

This way we make sure that when we implement actually another type of limiter, we will make sure that all methods are implemtend too.

@destogl sorry that I didn't leave any proper description in the PR. I went through the math inside your JointStaturationLimiter it is very well done for trajectories but the same cannot be applied to the CommandInterfaces and StateInterfaces

  • For instance, When you are in position control may be the velocity control is not active, then the desired velocity inside this handle will be zero and then basically you will make the position not move at all and also there are different cases that doesn't correspond to individual usecases. Likewise, there are other couple of things that mightn't work, so we will need one more thing for sure.
  • You are checking the dynamics constraints between the points, which is completely makes sense for those trajectories, and for the joint commands, we will have many issues. We can discuss about this.
  • We have to keep the joints data separate in the ResourceManager as if the joints belong to different HW components, the activation and deactivation of those particular joints shouldn't hinder the JointLimits in any way, so in this way it is more detached and modular in my opinion

What do you think about it?

@saikishor
Copy link
Author

@destogl thanks for taking time to do the review. I have left my comments, we can discuss it over here or over a call as you prefer.

@saikishor
Copy link
Author

saikishor commented Apr 15, 2024

After the call, We have decided to the merge the joint_range_limiter into the joint_saturation_limiter. So the idea is to reuse the header of the JointSaturationLimiter and create different .cpp files to have different plugin types, and this way we will be able to change the type and create plugins.

We have also discussed about adding the hard limits into the SoftLimits struct or create a whole new structure with hard_limits and optional soft limits, some thing like below

// We could think of a proper naming
struct JointURDFLimits
{
   std::optional<JointLimits> hard_limits_;
   std::optional<SoftJointLimits> soft_limits_;
}

@saikishor saikishor force-pushed the add/hw_joint_limiter branch from f1d5209 to cb115c6 Compare April 16, 2024 21:46
saikishor pushed a commit that referenced this pull request May 6, 2024
…r) (#6)

* Merge error handling possilibity on read and write.

* Ros2 control extensions rolling joint limits plugins (#5)

* Added initial structures for joint-limit plugins.

* Move Ruckig limiter to package joint_limits_enforcement_plugins and make it working.

Co-authored-by: AndyZe <zelenak@picknik.ai>

* Add option to automatically update parameters after getting them from parameter server.

* Modify simple joint limiting plugin (same as changes to moveit2 filter)

* Add backward_ros dependency for crash stack trace

* Check for required inputs in simple joint limiter

* Change services history QOS to 'keep all' so client req are not dropped

* Add missing on 'pluginlib' dependency explicitly.

* Update ControllerParameters structure to support custom prefix and use in filters.

* Update messge.

* Change controller param changed msg log level to info instead of error

---------

Co-authored-by: Denis Štogl <destogl@users.noreply.github.com>
Co-authored-by: AndyZe <zelenak@picknik.ai>
Co-authored-by: bijoua <bijou.abraham@technipfmc.com>
Co-authored-by: bijoua29 <73511637+bijoua29@users.noreply.github.com>
@saikishor saikishor force-pushed the add-simple-joint-limiter branch from 73dd1e1 to 3b3dcb3 Compare May 6, 2024 06:53
saikishor added 22 commits May 6, 2024 09:24
…uration limiter + merge them into a single library
@saikishor saikishor force-pushed the add/hw_joint_limiter branch from eee94bd to 415ea20 Compare May 6, 2024 07:28
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants